Skip to content

[Rough Locomotion] Part 2: H1/Cassie bipeds on Newton#5298

Open
hujc7 wants to merge 29 commits intoisaac-sim:developfrom
hujc7:jichuanh/rough-terrain-bipeds
Open

[Rough Locomotion] Part 2: H1/Cassie bipeds on Newton#5298
hujc7 wants to merge 29 commits intoisaac-sim:developfrom
hujc7:jichuanh/rough-terrain-bipeds

Conversation

@hujc7
Copy link
Copy Markdown

@hujc7 hujc7 commented Apr 16, 2026

1. Summary

Enable H1 and Cassie rough terrain on Newton by bumping the Newton pin,
upgrading mujoco-warp to 3.6.0, and restoring biped-specific reset
overrides that were lost in the parent PR's consolidation.

Chained on #5248 and #5289.

2. PhysX/Newton parity (1500 iter, 4096 envs, last30 avg)

Robot PhysX 1500 Newton 1500 Newton/PhysX
H1 +18.15 +24.05 132%
Cassie +19.57 +24.75 127%

Both bipeds in this PR reach parity or better on Newton at full 1500-iter
training. (300-iter smoke test results were misleading — Cassie read as 43%
at 300 iter but crossed PhysX decisively by 1500.)

3. h1 @ 3000-iter default (this PR ships h1's own max_iterations=3000)

The parity table above is from 1500-iter runs. h1's H1RoughPPORunnerCfg sets
max_iterations=3000 by default; re-running at that full iteration count confirms
and strengthens the Newton parity conclusion.

Backend r @ iter 2999 episode length ratio vs PhysX
Newton +26.83 1000.00 134%
PhysX +20.03 986.77 100%

Newton episode length pegged at 1000.00 (the env's episode_length_s upper bound)
= policy survives every full episode on every env — strong convergence signal.

3.1 Training curve (h1 on both backends)

iter Newton r / ep PhysX r / ep
300 11.29 / 983 7.86 / 922
500 13.68 / 957 4.00 / 938
1000 19.16 / 976 10.18 / 995
1500 24.54 / 993 16.98 / 982
2000 26.14 / 998 18.10 / 979
2500 26.83 / 1000 20.41 / 994
2999 26.83 / 1000 20.03 / 987

Newton reaches PhysX's iter-3000 final reward (20.03) by iter 1000 and plateaus
at 26.83 by iter 2500. PhysX is still climbing at iter 3000.

4. Newton pin bump: 2684d75381781c2 (1.1.0.dev0 → 1.2.0.dev0)

Needed. On pinned Newton 1.1.0, both bipeds in this PR fail regardless
of tuning (H1 = −5.75, Cassie = −4.62 at 300 iter). Bumping Newton enables
biped training; the exact commit responsible hasn't been bisected.

The range 2684d75..381781c2 spans 42 commits. Combined with the
default_shape_margin fix introduced in the parent chain (#5289 +
#5248's shared RoughPhysicsCfg), the bipeds now train. Both the margin
fix and the version bump contribute; attributing the win to either alone
is unverified.

Notable candidate commits in the bump range:

4.1 Breaking API changes in 1.2.0 (verified non-blocking)

All quadrupeds (Go1, Go2, A1, Anymal-B/C) and H1/Cassie pass on 1.2.0:

  • rigid_contact_normal standardized to A→B direction
  • body_qd realigned to COM-referenced linear velocity
  • shape_heightfield_datashape_heightfield_index / heightfield_data
  • SensorContact: include_totalmeasure_total
  • wp.array(dtype=X)wp.array[X] syntax

5. mujoco-warp dependency bump: 3.5.0.2 → 3.6.0

Newton 381781c2 depends on mujoco-warp~=3.6.0. Installing Newton with
--no-deps leaves an older mujoco-warp in place, causing
WarpCodegenKeyError: 'mjc_body_to_newton' undefined on biped init. The
setup.py in source/isaaclab_newton already pulls 3.6.0 transitively;
mentioning here because the --no-deps install path is a known foot-gun
during env maintenance.

6. Per-biped changes

Restore reset_robot_joints.params["position_range"] = (1.0, 1.0) for the
bipeds. Parent PR's event consolidation (07265de5f17) dropped these
overrides, causing the base default (0.5, 1.5) to scale precise biped init
poses by 50–150% on every reset — breaking the init state.

  • H1: restore position_range=(1.0, 1.0)
  • Cassie: restore position_range=(1.0, 1.0) + add
    actuators["legs"].armature=0.02 Newton-only preset for stability

7. Re-enable add_base_mass on H1 and Cassie

Both bipeds previously had self.events.add_base_mass = None — a pre-existing
convention from 2024-06 (PR #444 initial H1 locomotion) that was never revisited
even though the underlying reason is specific to each robot. With the parent
PR #5248 switching the shared default to log-uniform scale (1/1.25, 1.25)
(scale-invariant, geometric mean 1.0), the randomization is safer across robot
sizes — ±25% on H1's 15 kg torso is much gentler than the old (-5, 5) kg
absolute range.

7.1 H1: inherits shared default

No override needed. H1 torso ≈ 15 kg; ±25% scale range (11-19 kg) well within
the controller's robustness margin. H1 reward at iter 1499 (Newton):

  • add_base_mass = None (prior): +23.58
  • log-uniform scale (this PR): +24.02 (1.02× — essentially equal)

7.2 Cassie: (1.0, 1.25) heavier-bias override

Cassie's closed-loop Achilles rod coupling + hip PD tuning destabilize on
lighter-than-nominal pelvis mass (lower inertia → higher angular
acceleration per torque → overshoot → fall). Restricting the distribution
to [1.0, 1.25] log-uniform — never lighter, up to +25% heavier — preserves
most of the randomization benefit while avoiding the failure mode.

Ablation (Cassie, 1500-iter Newton, 4096 envs, seed 42):

Variant reward ep len vs None
None (prior default) 23.93 910 1.00×
(1/1.25, 1.25) sym25 14.15 850 0.59× ❌
(1/1.10, 1.10) tight10 14.53 831 0.61× ❌
(1.0, 1.25) heavier25 21.50 932 0.90×

Tightening the range symmetrically (tight10 ≈ sym25) did not help — the
magnitude isn't the issue, the lighter side is. Episode length actually
increases with randomization (932 vs 910 disabled), meaning the policy
is more stable during episodes — the lower aggregate reward is the
regularizer tax (more dof_torques_l2 paid handling heavier instances),
not degraded task completion.

8. Out of scope (separate follow-up PRs)

G1 and Digit are not in this PR's scope. Both require additional
tuning and/or upstream Newton work; moving them out of this PR so
H1/Cassie can merge independently.

  • G1 follow-up → tracked as WIP in [WIP][Rough Locomotion] Part 3: G1 on Newton (max_iterations 3000→5000, no physics tuning) #5312. Summary of findings:
    Removing 14 finger joints from the action space takes G1 PhysX from
    +11.68 → +20.54 (trains cleanly, beats H1 PhysX). G1 Newton still lags
    at ~47% of PhysX after Newton-only armature + damping presets; residual
    gap is physics-level and needs deeper work.
  • Digit: reward-shape overpenalization on PhysX is tractable (disabling
    lin_vel_z_l2 + removing stand_still / no_jumps lifts +0.80 → +14.22)
    but out of scope here. Digit Newton has a structural issue — digit_v4.usd
    contains connect equality constraints but they don't appear to be loaded
    by Newton's USD → Model importer, leaving 38 closed-loop DoFs free.
    Robot falls within 9 sim steps on every episode. Tracking separately; no
    config knob closes this gap.

The position_range=(1.0, 1.0) restore is still applied to G1 and Digit in
this PR as a minimal init-state sanity fix (the base-default scaling is an
unambiguous regression from parent PR #5248), but no training-quality claim
is made for those robots here.

9. Test plan

  • H1 300-iter Newton 1.2.0: reward +12.78 (beats PhysX +6.89) ✓
  • H1 1500-iter Newton 1.2.0: reward +24.05, 132% of PhysX ✓
  • Cassie 300-iter Newton 1.2.0: reward +6.11 (undersells 1500-iter ceiling)
  • Cassie 1500-iter Newton 1.2.0: reward +24.75, 127% of PhysX ✓
  • All quadruped results from [Rough Locomotion] Part 1: Quadrupeds on Newton #5248 unchanged on 1.2.0

10. Dependencies

ooctipus and others added 23 commits April 9, 2026 14:00
The ShapeConfig field is ``margin``, not ``contact_margin``. The
incorrect name silently created a dead attribute so the intended 1 cm
default shape margin was never applied, degrading contact quality on
triangle-mesh terrain for lightweight robots.
Consolidate per-env Newton solver settings into a shared RoughPhysicsCfg
in the base LocomotionVelocityRoughEnvCfg, removing duplicated config
from each robot's rough_env_cfg.

Per-robot overrides:
- Go1: armature=0.02 Newton preset for training stability
- Go2: njmax=400/nconmax=200 to prevent constraint budget overflow
- All non-"base" robots: body name overrides for base_com event

Also adds a Hydra preset regression test for the Go1 armature config.
@github-actions github-actions Bot added the documentation Improvements or additions to documentation label Apr 16, 2026
@github-actions github-actions Bot added the isaac-mimic Related to Isaac Mimic team label Apr 16, 2026
@greptile-apps
Copy link
Copy Markdown
Contributor

greptile-apps Bot commented Apr 16, 2026

Greptile Summary

This PR enables H1 and Cassie rough-terrain training on Newton by bumping the Newton pin to 1.2.0.dev0, restoring biped position_range=(1.0,1.0) resets lost in the parent consolidation, re-enabling add_base_mass randomization with an asymmetric (1.0,1.25) distribution for Cassie, and refactoring all robot configs to use inline __post_init__ overrides instead of the PresetCfg subclass pattern.

  • P1 — install conflict: setup.py pins mujoco-warp==3.5.0.2 while Newton 1.2.0.dev0 requires mujoco-warp~=3.6.0; pip's modern resolver will raise ResolutionImpossible on pip install -e \".[all]\".
  • P1 — runtime crash on PhysX: body_lin_vel_out_of_limit (and body_ang_vel_out_of_limit) call wp.to_torch() on asset.data.body_lin_vel_w, which is already a torch.Tensor on the PhysX backend — wp.to_torch() only accepts Warp arrays and will raise TypeError on every PhysX training run.

Confidence Score: 3/5

Not safe to merge: two P1 defects (mujoco-warp version conflict breaking installation, and wp.to_torch misuse crashing PhysX runs) must be resolved first.

Two independent P1 issues: the mujoco-warp pin conflict makes the newton extras uninstallable via standard pip, and the wp.to_torch() call in the core terminations file crashes every PhysX-backend training run that reaches the body velocity termination check. Both are on the changed code path with clear failure conditions.

source/isaaclab_newton/setup.py (mujoco-warp version conflict) and source/isaaclab/isaaclab/envs/mdp/terminations.py (wp.to_torch on torch tensor)

Important Files Changed

Filename Overview
source/isaaclab_newton/setup.py Newton pin bumped to 381781c2 (1.2.0.dev0) but mujoco-warp is still pinned to 3.5.0.2, conflicting with Newton 1.2.0's ~=3.6.0 requirement; also uses abbreviated commit SHA.
source/isaaclab/isaaclab/envs/mdp/terminations.py Adds body_lin_vel_out_of_limit and body_ang_vel_out_of_limit using wp.to_torch() on asset data that is a plain torch.Tensor on PhysX — will raise TypeError on every PhysX run.
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py Consolidates startup events into base EventsCfg, introduces shared RoughPhysicsCfg, adds body_lin_vel termination, and sets default events=EventsCfg() in LocomotionVelocityRoughEnvCfg.
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/h1/rough_env_cfg.py Restores position_range=(1.0,1.0) and correct base-body overrides for H1; removes old PresetCfg pattern in favor of inline post_init configuration.
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/cassie/rough_env_cfg.py Restores position_range=(1.0,1.0), adds Newton-only armature preset, sets asymmetric (1.0,1.25) mass randomization; stray double blank line.
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py Removes PresetCfg pattern; restores position_range=(1.0,1.0) and correct base-body event overrides for G1.
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py Removes PresetCfg pattern; adds explicit actuator joint list to fix 74 vs 64 DoF mismatch; out-of-scope for Newton parity claim.
source/isaaclab_newton/docs/CHANGELOG.rst Adds 0.5.15 entry documenting the Newton pin bump and mujoco-warp 3.6.0 dependency; version jumps from 0.5.13 to 0.5.15 matching extension.toml.

Flowchart

%%{init: {'theme': 'neutral'}}%%
flowchart TD
    A[LocomotionVelocityRoughEnvCfg] -->|inherits| B[EventsCfg\n physics_material\n add_base_mass body=base\n base_com preset newton=None\n collider_offsets\n reset_robot_joints]
    A -->|sim| C[RoughPhysicsCfg\n PhysX: gpu_max_rigid_patch_count\n Newton: MJWarpSolverCfg]

    B --> D[H1RoughEnvCfg\n body=torso_link\n position_range=1,1\n base_com=None]
    B --> E[CassieRoughEnvCfg\n body=pelvis\n position_range=1,1\n mass 1.0-1.25\n armature preset newton=0.02]
    B --> F[G1RoughEnvCfg\n body=torso_link\n add_base_mass=None\n position_range=1,1]
    B --> G[Go1/Go2RoughEnvCfg\n body=trunk/base\n armature preset newton=0.02]
    B --> H[A1/AnymalB/C/D\n body override per robot]

    A --> I[TerminationsCfg\n body_lin_vel_out_of_limit\n max_velocity=20 m/s]
    I -->|wp.to_torch P1| J{{Crash on PhysX:\nbody_lin_vel_w is\nalready torch.Tensor}}
Loading

Reviews (2): Last reviewed commit: "Re-enable add_base_mass on H1/Cassie wit..." | Re-trigger Greptile

# scene
self.scene.robot = CASSIE_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# Cassie armature for biped stability on rough terrain
self.scene.robot.actuators["legs"].armature = 0.02
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

P1 Armature applied to all backends, not Newton-only

actuators["legs"].armature = 0.02 is set unconditionally, so it also modifies the PhysX backend's Cassie env. Every other robot that uses a backend-specific armature (Go1, AnymalC) wraps the value in preset(default=0.0, newton=0.02, physx=0.0). If this is intentional for PhysX too, a comment explaining why would help; if it's Newton-only, it should use a preset to avoid silently changing the existing PhysX training baseline.

Suggested change
self.scene.robot.actuators["legs"].armature = 0.02
self.scene.robot.actuators["legs"].armature = preset(default=0.0, newton=0.02, physx=0.0)

^^^^^

* Added Newton rough terrain support for all remaining locomotion velocity
envs (Go1, Go2, A1, H1, Cassie, Anymal-B/C, G1, Digit).
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

P1 CHANGELOG overstates G1/Digit Newton support

The entry says Newton rough terrain is added for G1 and Digit, but the PR description documents that both still fail on the current Newton build (G1: ep_len=899 / reward=-6.97; Digit: ep_len=7 / reward=-3.25) due to pre-existing config issues. Including them in an "Added" bullet misleads users into thinking those envs are ready. Consider revising the bullet to only credit H1 and Cassie, and add a note for G1/Digit as a known issue.

Comment on lines 1 to +14
Changelog
---------

0.5.14 (2026-04-16)
~~~~~~~~~~~~~~~~~~~

Fixed
^^^^^

* Fixed incorrect attribute name ``contact_margin`` on Newton
``ShapeConfig`` in
:meth:`~isaaclab_newton.physics.NewtonManager.create_builder`. The
correct field is ``margin``. The typo created a dead attribute so the
intended 1 cm default shape margin was never applied.
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

P2 Missing CHANGELOG entry for Newton pin bump

setup.py bumps the Newton dependency from commit 2684d75 (1.1.0.dev0) to 381781c2 (1.2.0.dev0), but the current isaaclab_newton changelog top entry (0.5.14) only documents the contact_margin typo fix. Per the project's guidelines, every source-directory change requires a new version heading and entry. The pin bump — particularly the breaking API changes it carries (rigid_contact_normal direction flip, body_qd realignment, shape_heightfield_data rename, SensorContact.measure_total, new wp.array[X] syntax) — warrants its own Changed section in a new 0.5.15 release.

hujc7 pushed a commit to hujc7/IsaacLab that referenced this pull request Apr 18, 2026
- Drop Go2 njmax/nconmax override claim (not in rough_env_cfg code).
- Narrow scope to quadrupeds; biped support is in follow-up PR isaac-sim#5298.
hujc7 added 2 commits April 18, 2026 10:27
- Drop Go2 njmax/nconmax override claim (not in rough_env_cfg code).
- Narrow scope to quadrupeds; biped support is in follow-up PR isaac-sim#5298.
Go2 Newton was training to +6.86 on 1500 iter vs +13.73 PhysX (50% parity).
Missing armature preset caused under-damped joint oscillation: dof_acc_l2 penalty
was -0.35 (vs Go1 -0.12), 30% base_contact terminations, terrain curriculum
stuck at 1.22.

Mirroring Go1's existing preset (armature=0.02 for newton, default 0.0) lifts
Go2 Newton to +18.58 on 1500 iter — 135% of PhysX baseline, 98% of Go1 Newton.
PhysX path unchanged.

Also drops the redundant 'physx=0.0' key from Go1's preset since it restates
the default. The preset is now Newton-only, consistent with convention.
Copy link
Copy Markdown

@isaaclab-review-bot isaaclab-review-bot Bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Code Review: PR #5298 — Enable H1/Cassie rough terrain on Newton (pin bump)

Thank you for this substantial PR that enables H1 and Cassie bipeds on rough terrain for Newton with an impressive +127-132% PhysX parity score! The new FrameView architecture is well-designed. Below is a detailed review covering correctness, simplicity, and completeness.


✅ What Looks Good

  1. FrameView Architecture — Clean abstract base class (BaseFrameView) with well-defined contracts and backend-specific implementations (USD, Fabric, Newton). The factory pattern in FrameView automatically selects the correct backend at runtime.

  2. Comprehensive Contract Tests — The test_frame_view_contract.py defines invariants that all backends must satisfy, with separate test files for each backend. This is excellent for ensuring parity.

  3. Newton GPU Kernels — The Warp kernels in NewtonSiteFrameView are correctly designed for GPU-resident pose computation with proper handling of world-attached sites (site_body == -1).

  4. Sensor Refactoring — The _resolve_and_spawn helper in sensor_base.py elegantly handles the physics-body-to-child-prim redirection with a clear behavior matrix documented in the docstring.

  5. New Terminations — The body_lin_vel_out_of_limit and body_ang_vel_out_of_limit terminations correctly check for NaN velocities (solver singularities) in addition to magnitude limits.

  6. Config Consolidation — Moving startup events into the base EventsCfg reduces duplication across robot configs and makes the preset system more maintainable.


🔶 Suggestions / Minor Issues

1. Deprecation Warning Removal for attach_yaw_only

The deprecation warning code for attach_yaw_only was removed from ray_caster.py, but the attribute definition and its docstring remain in ray_caster_cfg.py. This leaves a deprecated attribute that now silently does nothing.

Suggestion: Either:

  • Keep the deprecation warning code to give users a migration path, OR
  • Remove the attribute entirely from RayCasterCfg (breaking change, but cleaner)
# In ray_caster_cfg.py — attribute still exists but is now a no-op:
attach_yaw_only: bool | None = None

2. Cassie-Specific Armature Setting

The armature adjustment for Cassie is applied directly to the actuator config:

# cassie/rough_env_cfg.py
self.scene.robot.actuators["legs"].armature = 0.02

This modifies the shared CASSIE_CFG object, which could leak to other configs if they reuse the same config instance.

Suggestion: Use .replace() or ensure CASSIE_CFG is always copied:

self.scene.robot = CASSIE_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# Then modify the copy

3. Test Coverage for _resolve_and_spawn

The new _resolve_and_spawn method in sensor_base.py has a well-documented behavior matrix, but I didn't see dedicated unit tests for all the documented paths (physics body redirect, non-physics existing prim, spawn at non-existing path, etc.).

Suggestion: Add unit tests covering each row of the behavior matrix to prevent regressions.

4. Potential Race Condition in FabricFrameView

In FabricFrameView.__init__, there's a physics event callback registration:

self._physics_event_callback = sim_ctx.physics_manager.subscribe_physics_event(...)

If the view is created after physics stepping has already begun, ensure the initial state is properly synchronized.


🔍 Questions for Clarification

  1. Breaking API Change: The removal of ray_cast_utils.py and _obtain_trackable_prim_view removes the automatic ArticulationView/RigidBodyView creation logic. Is this intentional? Users who relied on this auto-detection will now need to update their code.

  2. Newton Collision Pipeline: The new NewtonCollisionPipelineCfg(max_triangle_pairs=2_500_000) is a significant memory allocation. Is this value empirically tuned for rough terrain, or should it be documented as a tuning parameter?

  3. PhysX Parity at Higher Iterations: The parity results show Newton at 127-132% of PhysX reward. Was this with matched solver iteration counts? It would be helpful to note if Newton required different solver settings to achieve stability.


📋 Checklist

  • Newton pin bump version verified (381781c2 → 1.2.0.dev0)
  • mujoco-warp version updated to 3.6.0
  • FrameView contract tests pass for all backends
  • Biped reset position_range fixed to (1.0, 1.0)
  • Documentation updated for new terminations
  • CI labeler check passes

Summary

This is a well-structured PR that successfully enables biped locomotion on rough terrain for Newton. The FrameView abstraction is a solid architectural improvement. The main suggestions are around cleaning up the deprecated attach_yaw_only attribute and adding test coverage for the new _resolve_and_spawn helper.

Recommendation: Approve with minor suggestions addressed.

The feet_slide change in 07265de added `asset_cfg.body_ids[:contacts.shape[1]]`
to work around an assumed Newton body-name duplication for closed-loop bodies.
Verified empirically: USD has 2 bodies matching `.*_leg_toe_roll` on both
backends; the regex does not over-match `.*_rod_roll` auxiliary joints. The
slicing was unnecessary and crashed with the default `SceneEntityCfg('robot')`
(where body_ids is `slice(None)`) — flagged by review bot.

Fixes:
- rewards.py: restore `body_lin_vel_w[:, asset_cfg.body_ids, :2]`
- digit/rough_env_cfg.py: restore regex `body_names='.*_leg_toe_roll'`
  matching the sensor_cfg pattern; remove misleading comment.

Tested: Digit PhysX 10-iter and Digit Newton 5-iter both run feet_slide
without crashes.
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-bipeds branch from 43520bc to 7f8a773 Compare April 20, 2026 10:24
@kellyguo11 kellyguo11 moved this to In review in Isaac Lab Apr 20, 2026
hujc7 added a commit to hujc7/IsaacLab that referenced this pull request Apr 22, 2026
…verrides)

Change EventsCfg.add_base_mass from additive (-5, 5) kg uniform to
multiplicative (1/1.25, 1.25) log-uniform scale with distribution="log_uniform"
and operation="scale". The range is symmetric in log space (geometric mean
= 1.0), so the randomization has no net mass bias and is scale-invariant
across robot sizes — a single default works for the 2 kg pelvis of Cassie
and the 32 kg base of Anymal-D without per-robot tuning.

Drop the per-robot (-1.0, 3.0) additive overrides on A1, Go1, Go2 (introduced
in PR isaac-sim#3308 [Newton] Locomotion Velocity-Flat envs, 2025-09-18) which have
a +1 kg mean shift that biases controllers toward always-heavier nominal —
a 10% bias on A1's 10 kg base that was actively hurting convergence.

## Why the change

The old (-5, 5) kg additive default was a reasonable tune for Anymal-D
(≈16% range) but too wide for A1 (≈50%) and too narrow for H1 (≈10%).
PR isaac-sim#3308 addressed this with per-robot (-1, 3) overrides on small quadrupeds,
but the range remained asymmetric (mean shifted +1 kg) and tuning was
per-robot.

A multiplicative scale is more physically meaningful — mass scales in
ratio with actuator torque and gravity response, so the perturbation's
effect on gait is a fixed fraction regardless of robot mass. Log-uniform
over [1/1.25, 1.25] gives symmetric perturbation in log space with
geometric mean = 1.0, so the training distribution is unbiased.

## Ablation results (1500-iter Newton unless noted)

| Robot       | old default | new log-uniform | Δ           |
|-------------|------------:|----------------:|------------:|
| A1 @300     |        3.25 |           10.00 |       3.08x |
| Go1 @300    |       16.30 |           22.29 |       1.37x |
| Anymal-B @300 |      10.92 |           12.47 |       1.14x |
| Anymal-C @300 |      12.31 |           14.64 |       1.19x |
| Go2 @1499   |       18.58 |           24.71 |       1.33x |
| Anymal-D @1499 |     15.62 |           16.09 |       1.03x |

A1's 3x gain is the bias-removal effect: the old (-1, 3) applied +10%
mean mass shift on a 10 kg robot, forcing the controller to spend capacity
compensating for a nonphysical average instead of learning the nominal
gait. The new default's geometric mean 1.0 removes that bias entirely.

Biped configurations (H1, Cassie) are handled in the follow-up PR isaac-sim#5298.
Cassie specifically requires an asymmetric heavier-bias override due to
its closed-loop Achilles coupling being mass-sensitive; that override
ships alongside the biped changes.
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-bipeds branch from 7f8a773 to 09e0418 Compare April 22, 2026 08:00
…verrides)

Change EventsCfg.add_base_mass from additive (-5, 5) kg uniform to
multiplicative (1/1.25, 1.25) log-uniform scale with distribution="log_uniform"
and operation="scale". The range is symmetric in log space (geometric mean
= 1.0), so the randomization has no net mass bias and is scale-invariant
across robot sizes — a single default works for the 2 kg pelvis of Cassie
and the 32 kg base of Anymal-D without per-robot tuning.

Drop the per-robot (-1.0, 3.0) additive overrides on A1, Go1, Go2 (introduced
in PR isaac-sim#3308 [Newton] Locomotion Velocity-Flat envs, 2025-09-18) which have
a +1 kg mean shift that biases controllers toward always-heavier nominal —
a 10% bias on A1's 10 kg base that was actively hurting convergence.

## Why the change

The old (-5, 5) kg additive default was a reasonable tune for Anymal-D
(≈16% range) but too wide for A1 (≈50%) and too narrow for H1 (≈10%).
PR isaac-sim#3308 addressed this with per-robot (-1, 3) overrides on small quadrupeds,
but the range remained asymmetric (mean shifted +1 kg) and tuning was
per-robot.

A multiplicative scale is more physically meaningful — mass scales in
ratio with actuator torque and gravity response, so the perturbation's
effect on gait is a fixed fraction regardless of robot mass. Log-uniform
over [1/1.25, 1.25] gives symmetric perturbation in log space with
geometric mean = 1.0, so the training distribution is unbiased.

## Ablation results (1500-iter Newton unless noted)

| Robot       | old default | new log-uniform | Δ           |
|-------------|------------:|----------------:|------------:|
| A1 @300     |        3.25 |           10.00 |       3.08x |
| Go1 @300    |       16.30 |           22.29 |       1.37x |
| Anymal-B @300 |      10.92 |           12.47 |       1.14x |
| Anymal-C @300 |      12.31 |           14.64 |       1.19x |
| Go2 @1499   |       18.58 |           24.71 |       1.33x |
| Anymal-D @1499 |     15.62 |           16.09 |       1.03x |

A1's 3x gain is the bias-removal effect: the old (-1, 3) applied +10%
mean mass shift on a 10 kg robot, forcing the controller to spend capacity
compensating for a nonphysical average instead of learning the nominal
gait. The new default's geometric mean 1.0 removes that bias entirely.

Biped configurations (H1, Cassie) are handled in the follow-up PR isaac-sim#5298.
Cassie specifically requires an asymmetric heavier-bias override due to
its closed-loop Achilles coupling being mass-sensitive; that override
ships alongside the biped changes.
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-bipeds branch from 09e0418 to bf724d2 Compare April 22, 2026 08:03
hujc7 added 2 commits April 22, 2026 08:03
Bump Newton pin from 2684d75 (1.1.0) to 381781c2 (1.2.0) to fix biped
contact quality on triangle-mesh terrain. H1 and Cassie fail on 1.1.0
but train on 1.2.0.

Per-biped fixes (restore overrides dropped in parent PR's consolidation):
- All bipeds (H1, Cassie, G1, Digit): restore
  reset_robot_joints.params["position_range"] = (1.0, 1.0) — bipeds have
  precise init poses that should not be randomly scaled.
- Cassie: add leg armature=0.02 for stability on rough terrain.

Out of scope (pre-existing config issues, fail on PhysX too):
- G1: barely trains on PhysX (reward=0.14, 300 iter) — finger joints
  in action space dilute learning. Needs separate PR.
- Digit: falls in 7 steps on both Newton and PhysX — closed-loop
  kinematics / init pose issue. Needs separate PR.
Restore base-mass randomization on H1 and Cassie that was disabled with
add_base_mass = None in their rough-terrain configs (pre-existing biped
convention from 2024-06 PR isaac-sim#444, later reinforced by PR isaac-sim#4165's Newton NaN
TODO). The parent PR isaac-sim#5248 switches the shared default to log-uniform scale
(1/1.25, 1.25), which is safer for bipeds than the old additive (-5, 5) kg
(effectively ±25% on H1's torso vs ±100% on Cassie's pelvis).

- H1 inherits the shared default (symmetric ±25% scale, body_names="torso_link").
- Cassie overrides to (1.0, 1.25) asymmetric heavier-bias: lighter-than-
  nominal pelvis destabilizes Cassie's closed-loop Achilles rod coupling
  and hip PD response, while heavier-than-nominal dampens dynamics.

| Variant                        | reward | ep len | vs disabled |
|--------------------------------|-------:|-------:|------------:|
| None (disabled, prior default) |  23.93 |    910 |     1.00x   |
| (1/1.25, 1.25) sym25           |  14.15 |    850 |     0.59x x |
| (1/1.10, 1.10) tight10         |  14.53 |    831 |     0.61x x |
| **(1.0, 1.25) heavier25**      | **21.50** | **932** | **0.90x** |

Tightening the range symmetrically did not help (tight10 ~ sym25) — the
lighter side is what destabilizes, not the magnitude. Restricting to
[1.0, 1.25] (never lighter, up to +25% heavier) preserves most of the
randomization benefit while avoiding the failure mode. Episode length
also improves (932 vs 910), indicating the randomized policy is actively
more stable during episodes — the lower aggregate reward comes from extra
dof-torque regularizer paid to handle heavier instances, not degraded
task completion.

H1's larger base mass (≈15 kg torso) means ±25% on the default scale
(11-19 kg range) is well within the controller's robustness margin. H1
reward at iter 1499: 24.02 with mass rand on vs 23.58 with it disabled
(1.02x, essentially equal). Re-enabling provides sim-to-real robustness
at negligible training cost.
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-bipeds branch from bf724d2 to a2998e5 Compare April 22, 2026 08:04
@hujc7
Copy link
Copy Markdown
Author

hujc7 commented Apr 22, 2026

@greptileai Review — please re-review the latest commits (log-uniform mass randomization on #5248; biped H1/Cassie re-enable on #5298). Thanks.

@hujc7 hujc7 changed the title Enable H1/Cassie rough terrain on Newton (pin bump) [Rough Locomotion] Part 2: H1/Cassie bipeds on Newton Apr 22, 2026
Comment on lines 46 to +48
"mujoco-warp==3.5.0.2",
"PyOpenGL-accelerate==3.1.10",
"newton @ git+https://github.com/newton-physics/newton.git@2684d75bfa4bb8b058a93b81c458a74b7701c997",
"newton @ git+https://github.com/newton-physics/newton.git@381781c2",
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

P1 mujoco-warp pin conflicts with Newton 1.2.0 requirement

setup.py still pins mujoco-warp==3.5.0.2 while Newton 381781c2 (1.2.0.dev0) declares mujoco-warp~=3.6.0 in its own pyproject.toml. pip's modern resolver will raise ResolutionImpossible when both constraints are active, causing pip install -e ".[all]" to fail outright. The --no-deps footgun the PR description mentions is a symptom of the same root conflict.

Suggested change
"mujoco-warp==3.5.0.2",
"PyOpenGL-accelerate==3.1.10",
"newton @ git+https://github.com/newton-physics/newton.git@2684d75bfa4bb8b058a93b81c458a74b7701c997",
"newton @ git+https://github.com/newton-physics/newton.git@381781c2",
"mujoco==3.5.0",
"mujoco-warp~=3.6.0",
"PyOpenGL-accelerate==3.1.10",
"newton @ git+https://github.com/newton-physics/newton.git@381781c2",

Comment on lines +161 to +162
asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
) -> torch.Tensor:
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

P1 wp.to_torch() breaks on PhysX where body_lin_vel_w is already a torch tensor

wp.to_torch() accepts only Warp arrays — it does not accept torch tensors. On the PhysX backend asset.data.body_lin_vel_w is a regular torch.Tensor, so wp.to_torch(tensor) raises a TypeError at runtime. The same pattern applies to body_ang_vel_out_of_limit below. Since this termination is wired into TerminationsCfg shared by all robots and all backends (velocity_env_cfg.py:body_lin_vel), every PhysX training run that hits this termination code path will crash.

Replace with a direct tensor slice:

    body_vel = asset.data.body_lin_vel_w[:, asset_cfg.body_ids]

Copy link
Copy Markdown

@isaaclab-review-bot isaaclab-review-bot Bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

🤖 Isaac Lab Review Bot

Summary

This PR enables H1 and Cassie bipeds on rough terrain with Newton backend (achieving 127-132% of PhysX reward at 1500 iterations), introduces the new FrameView architecture with backend-agnostic pose queries, and re-enables base-mass randomization on bipeds with appropriate overrides. The implementation is solid with comprehensive training parity data.

Architecture Impact

FrameView refactoring: The new FrameView factory pattern (BaseFrameViewUsdFrameView, FabricFrameView, NewtonSiteFrameView) is a significant architectural improvement. The XformPrimView alias maintains backward compatibility. Multiple callers updated: isaaclab_mimic, terrain tests, ray caster sensors, interactive scene.

Biped config changes: H1 and Cassie now inherit from the consolidated EventsCfg base with log-uniform mass randomization. The position_range=(1.0, 1.0) fix for biped init poses is applied to all four bipeds (H1, Cassie, G1, Digit).

Cross-module impact: Low risk — changes are additive (new terminations, new FrameView backends) or consolidating existing patterns (mass randomization). The Newton pin bump (1.1.0 → 1.2.0) is required but API-compatible per the CHANGELOG notes.

Implementation Verdict

Ship it with conflict resolution — Clean implementation with well-documented training results. The FrameView architecture is well-designed with proper contract tests. The biped-specific overrides (Cassie armature, asymmetric mass randomization) are backed by empirical ablation data.

Test Coverage

Contract tests: test_frame_view_contract.py defines invariants all backends must satisfy (world/local pose consistency, indexed operations, parent-child relationships). Each backend (USD, Fabric, Newton) has its own test file importing these shared tests.

New terminations: body_lin_vel_out_of_limit and body_ang_vel_out_of_limit correctly check for NaN velocities (solver singularities) in addition to magnitude limits.

Hydra preset test: The existing test_hydra.py now tests the Go1 armature Newton preset.

🟡 Missing: The new _resolve_and_spawn helper in sensor_base.py has a well-documented behavior matrix but no dedicated unit tests covering all paths (physics body redirect, non-physics existing prim, spawn at non-existing path).

CI Status

  • labeler: ✅ pass
  • pre-commit/Build and Test: Not shown — may be pending or running on a different workflow

Branch Status

⚠️ This branch has merge conflicts (CONFLICTING / DIRTY merge state). The PR cannot be merged until conflicts are resolved. The author should rebase or merge from develop to resolve.

Findings

🔵 Improvement: source/isaaclab/isaaclab/sensors/sensor_base.py — Missing test coverage for _resolve_and_spawn
The new helper has a 5-row behavior matrix documented in the docstring, but no dedicated unit tests. Consider adding tests for each documented path to prevent regressions.

🟢 Note: Cassie armature applied directly to CASSIE_CFG.actuators
In cassie/rough_env_cfg.py:

self.scene.robot.actuators["legs"].armature = preset(default=0.0, newton=0.02)

This modifies the actuator config on the replaced robot config. Since CASSIE_CFG.replace() returns a copy and preset() creates a new PresetCfg, this is safe. No action needed.

🟢 Note: G1 disables mass randomization entirely
G1 sets self.events.add_base_mass = None while H1 uses the shared default and Cassie uses an asymmetric override. This is appropriate per the PR description (G1 needs separate tuning work tracked in #5312).

🟢 Note: Digit base_com references .default attribute

self.events.base_com.default.params["asset_cfg"].body_names = "torso_base"

This works because base_com is a PresetCfg with default=EventTerm(...), newton=None. Accessing .default is intentional to modify the PhysX-only event. Correct.


Recommendation: Resolve merge conflicts and this is ready to ship. The previous review's suggestions (deprecation warning for attach_yaw_only, test coverage for _resolve_and_spawn) remain valid but are minor improvements, not blockers.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

documentation Improvements or additions to documentation isaac-mimic Related to Isaac Mimic team

Projects

Status: In review

Development

Successfully merging this pull request may close these issues.

3 participants